SLAM User Guide

1. Configuration

Configuration file lies in config/ directory, stored in yaml format. Before you run the code, make sure you have correctly set the parameters.

  • 1.1 Sensor
    • imu: set to 0 means ignores IMU input, 1 means uses IMU input.

    • ins: set to 0 means ignores INSPVA input, 1 means uses INSPVA input.

    • num_of_cam: set to 1 means uses monocular camera, 2 means uses stereo camera.

    • cubicle: set to 0 means ignores object detection input, 1 means uses object detection input.

      Warning

      cubicle = 1 requires Cubicle Detection package to run meanwhile.

    • gps_initial: set to 1, then the initial robot body pose is aligned with GPS pose at the initial moment, for visualization and evaluation; otherwise SLAM starts at local frame.

    • imu_topic: set IMU topic name if use IMU data. IMU message is: sensor_msgs/Imu.

    • ins_topic: set INS topic name if use INS data. INSPVA message is: msg_novatel_inspva.

    • image0_topic: set left image topic name.

    • image1_topic: set right image topic name, if use stereo camera.

    • cubicle_topic: set object detection topic name, if enable cubicle flag. Cubicle message is: obstacle_msgs/MapInfo.

    • gps_topic: set GPS pose topic name, if enable gps_initial flag. GPS message has format geometry_msgs/PoseWithCovarianceStamped.

  • 1.2 Camera Calibration
    • estimate_extrinsic: set extrinsic parameter between IMU/INS and camera.

    • body_T_cam0: set extrinsic matrix from left camera to IMU/INS.

    • body_T_cam1: set extrinsic matrix from right camera to IMU/INS.

  • 1.3 Feature Extraction
    • use_gpu: set to 0 means use CPU to extract features; set to 1 means use GPU to accelerate.

    • use_gpu_acc_flow: set to 0 means use CPU to calculate optical flow; set to 1 means use GPU to accelerate.

      Note

      The above two settings set to 1 requires OpenCV installation with CUDA support. If you use native ROS OpenCV, there will be errors.

    • max_cnt: max feature number in feature tracking.

    • min_dis: minimal distance between two features.

    • F_threshold: RANSAC threshold based on fundamental matrix estimation.

  • 1.4 SLAM System Setting
    • multiple_thread: set to 1 means use multiple threading. 0 mode might be useful for debugging.

    • show_track: set to 1 means publish SLAM feature tracking image as a ROS image topic.

    • flow_back: set to 1 to perform forward and backward optical flow to improve feature tracking accuracy; set to 0 to save more time during tracking.

    • estimated_td: online optimization for the time offset between camera and IMU/INS.

    • td: initial value of time offset. unit: second. reading image clock + td = real image clock (IMU clock)

  • 1.5 Map Save & Load
    • load_previous_pose_graph: set to 1 means load and reuse prvious pose graph.

    • pose_graph_save_name: the path and map name to save to or load from.

2. Launch File

ROS Launch file lies in launch/ directory.

Note

If you play a ROS bag, please make the value of use_sim_time as true; otherwise, if you run live, please change it to false.

3. Demo on bus

  • If you want to run SSLAM solely, without the support of dynamic object filtering

    change cubicle in config file to 0 and run:

    roslaunch sslam_estimator bus.launch
    
  • If you want to run SSLAM Localization and Cubicle Detection together

    change cubicle in config file to 1 and run:

    roslaunch cubicle_detect demo.launch
    
  • Save Map

    In the terminal that is running SSLAM, type s then enter, a new map will be saved in the output folder.

  • Terminate the program

    In the terminal that is running SSLAM, type ctrl and c at the same time, the program will be shut down and the trajectory called vio.txt (SLAM realtime output) and vio_loop.txt (SLAM + loop closure + prior map optimization) are saved in output folder, together with gps.txt. Then you can use them to evaluate performance.

    Tip

    In the terminal that is running SSLAM, type n then enter, you will reset the program, and a new sequence will display from the point you reset it.

4. Demo on bus with GPS fusion

  • If you want to run SSLAM solely, without the support of dynamic object filtering

    change cubicle in config file to 0 and run:

    roslaunch sslam_estimator bus_global.launch
    
  • If you want to run SSLAM Localization and Cubicle Detection together

    change cubicle in config file to 1; change from bus_core.launch to bus_global_core.launch. Run:

    roslaunch cubicle_detect demo.launch
    
  • Save Map

    Same as section 3.

  • Terminate the program

    Same as section 3.

5. Visualization on OpenStreetMap

Clone the package ROS_leaflet_gps to a folder other than your catkin workspace.

  • Code Structure
    ROS_leaflet_gps
            ├── index.html                  # HTML front page
            ├── launch
            │   ├── LICENSE
            │   ├── novatel_fix.launch
            │   ├── novatel_opt.launch
            │   ├── novatel_pose.launch
            │   └── novatel_reuse.launch    # launch file to run with SSLAM
            ├── lib                         # Leaflet JS library for displaying map content
            ├── README.md
            ├── script_fix.js
            ├── scripts_opt.js
            ├── scripts_pose.js
            ├── scripts_resuse.js
            └── scripts_resuse_path.js      # JS script for our use
    
  • Open ROS Bridge Websocket to make Leaflet subscribe ROS messages
    roslaunch novatel_reuse.launch
    
  • Open OpenStreetMap to visualize trajectories

    Use internet explorer to open ROS_leaflet_gps/index.html.

6. Evaluation of SLAM results

  • Files to evaluate

    To evaluate the SLAM performance, find the 'TUM' format trajectory files vio_loop.txt and gps.txt in /output/ folder.

  • Evaluation Tool

    Install the package evo and follow the Wiki of evo to

evaluate in 'TUM' format.

  • Examples 1 - Evaluate Absolute Pose Error (ape) of Translation (unit: meter)

    . code-block:: bash

    mkdir stats evo_ape tum gps.txt vio_loop.txt -va –plot –plot_mode xy –save_results stats/soon_lee_Jun6_trans.zip

  • Examples 2 - Evaluate Relative Pose Error (rpe) of Rotation (unit: degree)

    . code-block:: bash

    mkdir stats evo_rpe tum gps.txt vio_loop.txt –pose_relation angle_deg –delta 1 –delta_unit m –plot –plot_mode xy –save_results stats/soon_lee_rot.zip